Note: This tutorial assumes that you have completed the previous tutorials: Multiple Tasks.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Wait on Multiple Tasks

Description: This tutorial shows you how to wait for all or any of a set of tasks.

Tutorial Level: BEGINNER

Next Tutorial: Wait on Conditions

Handling multiple tasks

In teer, most functions exist in versions taking multiple a list of task identifiers as input. In general, these function iterator apply the single-task version to every element of the list. However, in the case of waiting on multiple tasks, this is not so simple: Indeed, there are various possible semantics for waiting on more than one task. Should we stop waiting when any task finishes, or when all tasks finish? Teer proposes these two options through yield WaitAnyTasks and yield WaitAllTasks.

Waiting for any task to finish

The following code shows an exemple of waiting for any task to finish. It is inspired by an example code in teer's distribution:

   1 #!/usr/bin/env python
   2 import roslib; roslib.load_manifest('teer_tutorials')
   3 import rospy
   4 from teer_ros import *
   5 
   6 def main_task():
   7     def printer(nr):
   8         counter = 0
   9         while counter < nr:
  10             sched.printd(str(counter) + ' (on ' + str(nr) + ')')
  11             yield WaitDuration(0.5)
  12             counter += 1
  13         sched.printd(str(sched.exit_waiting))
  14 
  15     id1 = sched.new_task(printer(5))
  16     id2 = sched.new_task(printer(10))
  17     ret = yield WaitAnyTasks([id1,id2])
  18     print ret
  19     sched.kill_tasks([id1,id2])
  20 
  21 rospy.init_node('teer_wait_multiple')
  22 sched = Scheduler()
  23 sched.new_task(main_task())
  24 sched.run()

In this code, the main task creates two printer tasks, one counting up to 5 and the other counting up to 10. A counting task ends when it has finished counting. Using WaitAnyTasks, the main tasks blocks until the first counting tasks finishes, and then kills the remaining task. Note that it is safe to kill an already-dead tasks.

Waiting for all tasks to finish

If in the above code we replace WaitAnyTasks by WaitAllTasks the main task will block until all tasks have finished counting.

Beside time and tasks, it is also possible to wait on conditions, as we will see in the next tutorial.

Wiki: executive_teer/Tutorials/Wait Multiple (last edited 2012-02-24 15:21:35 by StephaneMagnenat)